-
Notifications
You must be signed in to change notification settings - Fork 91
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
[WIP] Testing of migration to ROS2 Humble #737
base: master
Are you sure you want to change the base?
Conversation
[558] FAILED on noeticdocker build failed |
template <typename T> | ||
void declare_dynamic_parameter(const std::string& name, T* const param, const T& default_value) |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
declare_dynamic_parameter()
function is added to replace dynamic_reconfigure
.
// This function is copied from the "jazzy" branch of rclcpp/src/rclcpp/node_interfaces/node_logging.cpp | ||
void NeonavigationNode::create_logger_services() |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
class TestTerminatingProcessStops(unittest.TestCase): | ||
|
||
def test_proc_terminates(self, proc_info: ActiveProcInfoHandler, test_cmd: Node) -> None: | ||
proc_info.assertWaitForShutdown( # type: ignore[no-untyped-call] | ||
process=test_cmd, timeout=120.0 | ||
) | ||
self.assertEqual(proc_info[test_cmd].returncode, 0) |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
This replaces the rostest. When test_safety_limiter
fails, it returns a value other than 0. This function waits for the test_safety_limiter
to finish and then checks the value returned.
set(ament_cmake_uncrustify_FOUND TRUE) | ||
set(ament_cmake_cpplint_FOUND TRUE) |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Currently, we are using clang-format, so these checks are disabled.
[559] FAILED on noeticdocker build failed |
, tfl_(tfbuf_) | ||
, last_cloud_stamp_(0, 0, get_clock()->get_clock_type()) |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
We need to use rclcpp::Time
carefully. It has a member variable named clock_type
, and comparing instances with different clock_types
throws an exception.
When an instance of the rclcpp::Time
class is contracted using the default constructor, clock_type
is RCL_SYSTEM_TIME. On the other hand, the clock_type of instances created by rclcpp::Node::now()
or by converting built_in_interfaces::msg::Time
is RCL_ROS_TIME.
Therefore, the following code throws an exception.
if (this->now() > rclcpp::Time())
To prevent this, it is necessary to explicitly set clock_type
in the constructor.
if (this->now() > rclcpp::Time(0, 0, get_clock()->get_clock_type()))
transform *= odom_to_path; | ||
transform_delay = (ros::Time::now() - transform.stamp_).toSec(); | ||
transform_delay = tf2::durationToSec(tf2_ros::fromRclcpp(now()) - transform.stamp_); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
In ROS2, the type of stamp_
of tf2::Stamped
is changed to tf2::TimePoint
. The conversion from tf2::TimePoint
to rclcpp::Time
should also be carefully performed.
The clock_type of the instance of rclcpp::Time
class created by tf2_ros::toRclcpp()
is RCL_SYSTEM_TIME, and an exception is thrown when compared to the instance created by rclcpp::Node::now()
.
Here, this problem is avoided by converting the return value of rclcpp::Node::now()
to tf2::TimePoint
.
const rclcpp::Time pcl_stamp = pcl_conversions::fromPCL(cloud_accum_->header.stamp); | ||
const bool can_transform = tfbuf_.canTransform(base_frame_id_, cloud_accum_->header.frame_id, pcl_stamp); | ||
const rclcpp::Time stamp = can_transform ? pcl_stamp : rclcpp::Time(0); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Note that the clock_type
of the instance created by pcl_conversions::fromPCL()
is also RCL_SYSTEM_TIME. Here, the problem does not occur because pcl_stamp
is only used as arguments for tf2 methods in which clock_type
is ignored.
[560] FAILED on noeticdocker build failed |
using std::chrono::duration_cast; | ||
using std::chrono::nanoseconds; | ||
|
||
class RosRate : public rclcpp::RateBase |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
rclcpp::Rate
ignores use_sim_time
option, so I added a new rate class to use the ROS-time clock.
Only trajectory_tracker and safety_limiter is updated.